Skip to content

Joystick improvements#14275

Open
AndKe wants to merge 1 commit intomavlink:masterfrom
AndKe:joystick
Open

Joystick improvements#14275
AndKe wants to merge 1 commit intomavlink:masterfrom
AndKe:joystick

Conversation

@AndKe
Copy link
Copy Markdown
Contributor

@AndKe AndKe commented Apr 10, 2026

Description

This solves #14274
1: Allows joysticks with "one way" axis, like "L2, R2" or playstation and other controllers, throttle sliders. if the user is unable to generate "opposite" input during calibration, the option is to click "unable".
2: This does not affect the standard 1-4 axis calibration, which still requires perfect input.
3: in advanced settings, there is a checkbox
image

This checkbox enables "RC_OVERRIDE" packets for the AUX channels.
This way, any payload can monitor RC_CHANNELS, and see not only MANUAL_CONTROL on ch 1-4 , but also the AUX channels (which are otherwise not emitted in the telemetry, and not observable by payload/companion computer)

Also: it solves

Type of Change

  • Bug fix (non-breaking change that fixes an issue)
  • New feature (non-breaking change that adds functionality)
  • Breaking change (fix or feature that would cause existing functionality to change)
  • Documentation update
  • Refactoring (no functional changes)
  • CI/Build changes
  • Other

Testing

  • Tested locally
  • Added/updated unit tests
  • Tested with simulator (SITL)
  • Tested with hardware

Platforms Tested

  • Linux
  • Windows
  • macOS
  • Android
  • iOS

Flight Stacks Tested

  • PX4
  • ArduPilot

Screenshots

Checklist

  • [x ] I have read the Contribution Guidelines
  • [ x] I have read the Code of Conduct
  • [ hopefully] My code follows the project's coding standards
  • I have added tests that prove my fix/feature works
  • New and existing unit tests pass locally

Related Issues


By submitting this pull request, I confirm that my contribution is made under the terms of the project's dual license (Apache 2.0 and GPL v3).

Copilot AI review requested due to automatic review settings April 10, 2026 17:40
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds support for “one-way” joystick axes during calibration (e.g., triggers/sliders) and introduces an optional mode to emit AUX1–AUX6 via RC_CHANNELS_OVERRIDE so companion/payload systems can observe AUX channel values.

Changes:

  • Adds an “Unable” button during optional extension low-step calibration to allow one-sided axis calibration.
  • Updates joystick axis normalization to handle one-sided calibrations and adds PWM mapping for AUX override output.
  • Adds a new joystick setting/UI toggle to enable RC_CHANNELS_OVERRIDE for AUX1–AUX6 and implements the vehicle-side message send/release behavior.

Reviewed changes

Copilot reviewed 12 out of 12 changed files in this pull request and generated 4 comments.

Show a summary per file
File Description
test/Joystick/JoystickTest.cc Extends unit coverage for one-sided axis normalization in _adjustRange.
src/Vehicle/VehicleSetup/RemoteControlCalibrationController.h Adds QML-facing API for “Unable” button visibility/click handling and optional-step skipping.
src/Vehicle/VehicleSetup/RemoteControlCalibrationController.cc Implements optional-step skip logic and validation adjustments for one-sided extension channels.
src/Vehicle/VehicleSetup/RemoteControlCalibration.qml Adds “Unable” button to the calibration UI, shown only on optional extension low steps.
src/Vehicle/VehicleSetup/JoystickComponentSettings.qml Adds advanced setting checkbox to enable AUX RC_CHANNELS_OVERRIDE.
src/Vehicle/Vehicle.h Adds new vehicle API for sending joystick AUX RC override data and tracks override active state.
src/Vehicle/Vehicle.cc Implements RC_CHANNELS_OVERRIDE send/release logic for AUX channels.
src/Settings/JoystickSettings.h Adds useRcOverrideForAuxChannels setting Fact.
src/Settings/JoystickSettings.cc Registers the new joystick setting Fact.
src/Settings/Joystick.SettingsGroup.json Defines metadata for the new setting (label/default).
src/Joystick/Joystick.h Adds helper declaration for mapping joystick axis values to RC override PWM.
src/Joystick/Joystick.cc Adds one-sided axis handling in _adjustRange, PWM conversion helper, and vehicle callout for AUX override.

Comment thread src/Joystick/Joystick.cc
Comment on lines +860 to +871
uint16_t Joystick::_adjustRangeToRcOverridePwm(int value, const AxisCalibration_t &calibration, bool withDeadbands)
{
const float normalizedValue = _adjustRange(value, calibration, withDeadbands);
const bool oneSidedAxis = (calibration.center == calibration.min) || (calibration.center == calibration.max);

float pwmValue = 1500.0f + (std::clamp(normalizedValue, -1.0f, 1.0f) * 500.0f);
if (oneSidedAxis) {
pwmValue = 1000.0f + (std::clamp(normalizedValue, 0.0f, 1.0f) * 1000.0f);
}

return static_cast<uint16_t>(std::lround(std::clamp(pwmValue, 1000.0f, 2000.0f)));
}
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_adjustRangeToRcOverridePwm uses std::lround, but this translation unit doesn’t include <cmath>. Depending on indirect includes, this can fail to compile (or compile inconsistently across platforms/compilers). Add the proper standard header for std::lround.

Copilot uses AI. Check for mistakes.
Comment thread src/Joystick/Joystick.cc
Comment on lines +860 to +871
uint16_t Joystick::_adjustRangeToRcOverridePwm(int value, const AxisCalibration_t &calibration, bool withDeadbands)
{
const float normalizedValue = _adjustRange(value, calibration, withDeadbands);
const bool oneSidedAxis = (calibration.center == calibration.min) || (calibration.center == calibration.max);

float pwmValue = 1500.0f + (std::clamp(normalizedValue, -1.0f, 1.0f) * 500.0f);
if (oneSidedAxis) {
pwmValue = 1000.0f + (std::clamp(normalizedValue, 0.0f, 1.0f) * 1000.0f);
}

return static_cast<uint16_t>(std::lround(std::clamp(pwmValue, 1000.0f, 2000.0f)));
}
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new PWM mapping path (_adjustRangeToRcOverridePwm) is untested. There are existing unit tests for _adjustRange, so it would be good to add tests that verify the 1000–2000µs mapping for both normal (-1..1) and one-sided (0..1) axes, including reversed calibration.

Copilot uses AI. Check for mistakes.
Comment thread src/Vehicle/Vehicle.cc
Comment on lines +4198 to +4202
0,
0,
static_cast<uint16_t>(UINT16_MAX - 1),
static_cast<uint16_t>(UINT16_MAX - 1),
0,
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The RC_CHANNELS_OVERRIDE packing uses UINT16_MAX - 1 (65534) for some “unused” channels (chan9/chan10), while other unused channels use 0. 65534 is not a standard MAVLink sentinel and is also far outside the valid 1000–2000µs PWM range, so if interpreted as an override it could produce an invalid command. Please use the MAVLink-defined ignore/release sentinel values consistently for all non-overridden channels (and consider using named constants to avoid mistakes).

Copilot uses AI. Check for mistakes.
Comment thread src/Vehicle/Vehicle.cc
Comment on lines +4231 to +4232
channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(UINT16_MAX - 1),
channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(UINT16_MAX - 1),
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same concern in the active override message: when Aux5/Aux6 are disabled, the code sends UINT16_MAX - 1 for chan9/chan10. Please verify the correct MAVLink sentinel for “ignore/release” on these fields and use it consistently (avoid 65534 unless the spec explicitly defines it).

Suggested change
channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(UINT16_MAX - 1),
channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(UINT16_MAX - 1),
channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(0),
channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(0),

Copilot uses AI. Check for mistakes.
@codecov
Copy link
Copy Markdown

codecov bot commented Apr 10, 2026

Codecov Report

❌ Patch coverage is 4.82759% with 138 lines in your changes missing coverage. Please review.
⚠️ Please upload report for BASE (master@77a19a4). Learn more about missing BASE report.

Files with missing lines Patch % Lines
...VehicleSetup/RemoteControlCalibrationController.cc 0.00% 53 Missing ⚠️
src/Joystick/Joystick.cc 13.46% 41 Missing and 4 partials ⚠️
src/Vehicle/Vehicle.cc 0.00% 39 Missing ⚠️
src/Settings/JoystickSettings.cc 0.00% 0 Missing and 1 partial ⚠️

❌ Your patch check has failed because the patch coverage (4.82%) is below the target coverage (30.00%). You can increase the patch coverage or adjust the target coverage.

Additional details and impacted files

Impacted file tree graph

@@            Coverage Diff            @@
##             master   #14275   +/-   ##
=========================================
  Coverage          ?   25.47%           
=========================================
  Files             ?      752           
  Lines             ?    68021           
  Branches          ?    31542           
=========================================
  Hits              ?    17327           
  Misses            ?    38074           
  Partials          ?    12620           
Flag Coverage Δ
unittests 25.47% <4.82%> (?)

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
src/Joystick/Joystick.h 15.55% <ø> (ø)
src/Vehicle/Vehicle.h 35.18% <ø> (ø)
.../VehicleSetup/RemoteControlCalibrationController.h 0.00% <ø> (ø)
src/Settings/JoystickSettings.cc 16.00% <0.00%> (ø)
src/Vehicle/Vehicle.cc 22.46% <0.00%> (ø)
src/Joystick/Joystick.cc 8.20% <13.46%> (ø)
...VehicleSetup/RemoteControlCalibrationController.cc 0.00% <0.00%> (ø)

Continue to review full report in Codecov by Sentry.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 77a19a4...3991cc3. Read the comment docs.

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.
  • 📦 JS Bundle Analysis: Save yourself from yourself by tracking and limiting bundle sizes in JS merges.

@github-actions
Copy link
Copy Markdown
Contributor

Build Results

Platform Status

Platform Status Details
Linux Passed View
Windows Passed View
MacOS Passed View
Android Passed View

All builds passed.

Pre-commit

Check Status Details
pre-commit Failed (non-blocking) View

Pre-commit hooks: 4 passed, 36 failed, 7 skipped.

Test Results

linux-coverage: 78 passed, 0 skipped
linux-sanitizers: 78 passed, 0 skipped
Total: 156 passed, 0 skipped

Code Coverage

Coverage: 58.0%

No baseline available for comparison

Artifact Sizes

Artifact Size
QGroundControl 247.82 MB
QGroundControl-aarch64 177.25 MB
QGroundControl-installer-AMD64 134.84 MB
QGroundControl-installer-AMD64-ARM64 77.45 MB
QGroundControl-installer-ARM64 106.18 MB
QGroundControl-linux 338.32 MB
QGroundControl-mac 188.81 MB
QGroundControl-windows 188.84 MB
QGroundControl-x86_64 172.36 MB
No baseline available for comparison

Updated: 2026-04-10 18:34:38 UTC • Triggered by: MacOS

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants